(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Adding a new detector to the recognition infrastructure

Description: This tutorial shows how to add a new detector to the recognition infrastructure

Keywords: rein, object detection

Tutorial Level: BEGINNER

Introduction

This tutorial show the process of adding a new object detector to the recognition pipeline. Check the recognition infrastructure wiki page to learn about the architecture of the pipeline.

In this tutorial we assume that we add a new object detection algorithm called 'Awesome' to the pipeline. When adding a new detector, two classes must be created: one that contains the algorithm and does all the heavy-lifting and a ROS nodelet that acts as a thin wrapper around the algorithm.

Start by going to the rein package:

roscd rein

Adding the object detector

The algorithm source will go into include/rein/algorithms/detection (the header file) and src/algorithms (the cpp file).

File include/rein/algorithms/detection/awesome_detector.h:

   1 #ifndef AWESOME_H_
   2 #define AWESOME_H_
   3 
   4 #include "rein/algorithms/detection/detector.h"
   5 
   6 namespace rein {
   7 
   8 class AwesomeDetector : public Detector
   9 {
  10 public:
  11     AwesomeDetector(ModelStoragePtr model_storage) : Detector(model_storage) {};
  12 
  13     /**
  14     * \brief Run the object detector.
  15     */
  16     virtual void detect();
  17 
  18     /**
  19     * Each detector will have an unique name. This returns the detector name.
  20     * @return name of the detector
  21     */
  22     virtual std::string getName() { return "Awesome"; }
  23 
  24     /**
  25     * Loads pre-trained models for a list of objects.
  26     * @param models list of objects to load
  27     */
  28     virtual void loadModels(const std::vector<std::string>& models);
  29 };
  30 }
  31 #endif /* AWESOME_H_ */
  32 

File src/algorithms/awesome_detector.cpp:

   1 #include <rein/algorithms/detection/awesome_detector.h>
   2 
   3 namespace rein
   4 {
   5 
   6 void AwesomeDetector::detect()
   7 {
   8     // Using the image_, point_cloud_ and masks_ fields as input data
   9     // and implement the 'awesome' object detection algorithm here
  10 
  11     // for example, you could use a sliding-window technique to search for
  12     // object in the current image
  13     int skip = 8;
  14     for (int y=0;y<image_.rows;y+=skip) {
  15         for (int x=0;x<image_.cols;x+=skip) {
  16             // look for object at image(x,y)
  17 
  18             // Store the resulting detections in the detections_ field.
  19             if (/*object found*/) {
  20                 Detection crt_detection;
  21                 crt_detection.label = /*object name*/;
  22                 crt_detection.mask.roi.x = x;
  23                 crt_detection.mask.roi.y = y;
  24                 crt_detection.mask.roi.width = /*object width*/;
  25                 crt_detection.mask.roi.height = /*object height*/;
  26                 crt_detection.score = /* confidence score */;
  27                 crt_detection.detector = getName();
  28 
  29                 detections_.detections.push_back(crt_detection);
  30             }
  31         }
  32     }
  33 }
  34 
  35 
  36 void AwesomeDetector::loadModels(const std::vector<std::string>& models)
  37 {
  38     for (size_t i=0;i<models.size();++i) {
  39         std::string model_blob;
  40         model_storage_->loadModel(models[i],getName(),model_blob);
  41 
  42         // the model is now stored in model_blob in some serialized form
  43         // it's the detector's job to serialize/deserialize the model
  44     }
  45 }
  46 
  47 }

The AwesomeDetector::detect() is the 'main' method of your detector, where all the work is done. It is assumed that when this method is called by the framework, the image_, point_cloud_ and masks_ fields of the base class have already be set to the correct values and they can be used by the detection algorithm. After the algorithm has finished processing the image/point cloud it should store the results in the detections_ field of the base class.

Adding the nodelet wrapper

The nodelet source will go into include/rein/nodelets (the header file) and src/nodelets (the cpp file).

File include/rein/nodelets/detection/awesome_nodelet.h:

   1 #ifndef AWESOME_NODELET_H_
   2 #define AWESOME_NODELET_H_
   3 
   4 #include "rein/nodelets/detection/detector.h"
   5 
   6 namespace rein {
   7 
   8 class AwesomeNodelet : public DetectorNodelet
   9 {
  10 public:
  11     /**
  12      * Initializes the nodelet
  13      */
  14     virtual void childInit(ros::NodeHandle& nh);
  15 };
  16 
  17 }
  18 #endif /* AWESOME_NODELET_H_ */
  19 

File src/nodelets/awesome_nodelet.cpp:

   1 #include "rein/nodelets/detection/awesome_nodelet.h"
   2 #include "rein/algorithms/detection/awesome_detector.h"
   3 #include "rein/algorithms/model_database.h"
   4 
   5 #include <pluginlib/class_list_macros.h>
   6 
   7 namespace rein
   8 {
   9 
  10 void AwesomeNodelet::childInit(ros::NodeHandle& nh)
  11 {
  12     use_image_ = true;
  13     use_point_cloud_ = false;
  14     use_masks_ = false;
  15 
  16     std::string db_type;
  17     nh.param<std::string>("db_type", db_type, "postgresql");
  18     std::string connection_string;
  19     if (!nh.getParam("connection_string", connection_string)) {
  20         ROS_ERROR("Parameter 'connection_string' is missing");
  21     }
  22     // instantiate the detector
  23     ModelStoragePtr model_storage = boost::make_shared<ModelDatabase>(db_type, connection_string);
  24     detector_ = boost::make_shared<AwesomeDetector>(model_storage);
  25 }
  26 
  27 }
  28 
  29 /**
  30 * Pluginlib declaration. This is needed for the nodelet to be dynamically loaded/unloaded
  31 */
  32 typedef rein::AwesomeNodelet AwesomeNodelet;
  33 PLUGINLIB_DECLARE_CLASS (rein, AwesomeNodelet, AwesomeNodelet, nodelet::Nodelet);

The above AwesomeNodelet class has only one method, childInit() where nodelet initialization code is placed. In the example above, for the 'Awesome' nodelet we set the default values for the use_image_, use_point_cloud_ and use_masks_ parameters, instructing the nodelet to only subscribe to images. These are only default values and can be overwritten at runtime using ROS parameters.

Next, we initialize the detector_ field with the type of detector we are wrapping (in this case rein::AwesomeDetector). The AwesomeDetector's constructor requires a ModelStorage implementation and for that we use the ModelDatabase object which can persist models to a database.

For the nodelet to be dynamically loaded/unloaded a PLUGINLIB_DECLARE_CLASS() macro must be added as in the example above. The nodelet class must be also included in the nodelet manifest file (in this case rein/nodelet.xml):

   1     <class name="rein/AwesomeNodelet" type="AwesomeNodelet" base_class_type="nodelet::Nodelet">
   2         <description>
   3             AwesomeNodelet runs an awesome object detector.
   4         </description>
   5     </class>

Launching the nodelet

The nodelet can be launched in standalone mode (mostly for debugging purposes), from the command line:

rosrun nodelet nodelet standalone rein/AwesomeNodelet __name:=awesome awesome/image:=/narrow_stereo/left/image_rect

or from a launch file:

   1 <launch>
   2     <node pkg="nodelet" type="nodelet" name="awesome" args="standalone rein/AwesomeNodelet" output="screen">
   3         <remap from="awesome/image" to="/narrow_stereo/left/image_rect" />
   4         <rosparam>
   5             db_type: postgresql
   6             connection_string: "host=wgs36 dbname=recognition_models user=willow password=willow"
   7         </rosparam>
   8     </node>
   9 </launch>

When using the detector on the robot it would be loaded together with other nodelets as part of the same process, using a nodelet manager (see the nodelet page for more details):

   1 <launch>
   2     <node pkg="nodelet" type="nodelet" name="rec_pipeline_manager" args="manager" output="screen" />
   3 
   4     <node pkg="nodelet" type="nodelet" name="awesome" args="load rein/AwesomeNodelet rec_pipeline_manager" output="screen">
   5         <remap from="awesome/image" to="/narrow_stereo/left/image_rect" />
   6         <rosparam>
   7             db_type: postgresql
   8             connection_string: "host=wgs36 dbname=recognition_models user=willow password=willow"
   9         </rosparam>
  10     </node>
  11 </launch>

Wiki: recognition_pipeline/Tutorials/Adding a new object detector in the recognition infrastructure (last edited 2011-03-23 10:08:35 by KoenBuys)